My Project
Loading...
Searching...
No Matches
JAKAZuRobot.h
1
8#ifndef _JAKAAPI_H_
9#define _JAKAAPI_H_
10
11#include <stdio.h>
12#include <string>
13#include <stdint.h>
14#include "jkerr.h"
15#include "jktypes.h"
16
17#if defined(_WIN32) || defined(WIN32)
21#if __cpluscplus
22
23#ifdef DLLEXPORT_API
24#undef DLLEXPORT_API
25#endif // DLLEXPORT_API
26
27#ifdef DLLEXPORT_EXPORTS
28#define DLLEXPORT_API __declspec(dllexport)
29#else // DLLEXPORT_EXPORTS
30#define DLLEXPORT_API __declspec(dllimport)
31#endif // DLLEXPORT_EXPORTS
32
33#else // __cpluscplus
34
35#define DLLEXPORT_API
36
37#endif // __cpluscplus
38
39#elif defined(__linux__)
40
41#define DLLEXPORT_API __attribute__((visibility("default")))
42
43#else
44
45#define DLLEXPORT_API
46
47#endif // defined(_WIN32) || defined(WIN32)
48
49class DLLEXPORT_API JAKAZuRobot
50{
51public:
56
62 errno_t login_in(const char *ip);
63
68 errno_t login_out();
69
74 errno_t power_on();
75
80 errno_t power_off();
81
86 errno_t shut_down();
87
92 errno_t enable_robot();
93
98 errno_t disable_robot();
99
109 errno_t jog(int aj_num, MoveMode move_mode, CoordType coord_type, double vel_cmd, double pos_cmd);
110
115 errno_t jog_stop(int num);
116
125 errno_t joint_move(const JointValue *joint_pos, MoveMode move_mode, BOOL is_block, double speed);
126
138 errno_t joint_move(const JointValue *joint_pos, MoveMode move_mode, BOOL is_block, double speed, double acc, double tol, const OptionalCond *option_cond);
139
148 errno_t linear_move(const CartesianPose *end_pos, MoveMode move_mode, BOOL is_block, double speed);
149
163 errno_t linear_move(const CartesianPose *end_pos, MoveMode move_mode, BOOL is_block, double speed, double accel, double tol, const OptionalCond *option_cond, double ori_vel=3.14, double ori_acc=12.56);
164
183 errno_t circular_move(const CartesianPose *end_pos, const CartesianPose *mid_pos, MoveMode move_mode, BOOL is_block, double speed, double accel, double tol, const OptionalCond *option_cond, int circle_cnt = 0, int circle_mode = 0);
184
190 errno_t servo_move_enable(BOOL enable);
191
198 errno_t servo_j(const JointValue *joint_pos, MoveMode move_mode);
199
207 errno_t servo_j(const JointValue *joint_pos, MoveMode move_mode, unsigned int step_num);
208
215 errno_t servo_p(const CartesianPose *cartesian_pose, MoveMode move_mode);
216
224 errno_t servo_p(const CartesianPose *cartesian_pose, MoveMode move_mode, unsigned int step_num);
225
233 errno_t set_digital_output(IOType type, int index, BOOL value);
234
242 errno_t set_analog_output(IOType type, int index, float value);
243
251 errno_t get_digital_input(IOType type, int index, BOOL *result);
252
260 errno_t get_digital_output(IOType type, int index, BOOL *result);
261
269 errno_t get_analog_input(IOType type, int index, float *result);
270
278 errno_t get_analog_output(IOType type, int index, float *result);
279
285 errno_t is_extio_running(BOOL *is_running);
286
291 errno_t program_run();
292
297 errno_t program_pause();
298
303 errno_t program_resume();
304
309 errno_t program_abort();
310
316 errno_t program_load(const char *file);
317
323 errno_t get_loaded_program(char *file);
324
330 errno_t get_current_line(int *curr_line);
331
337 errno_t get_program_state(ProgramState *status);
338
344 errno_t set_rapidrate(double rapid_rate);
345
351 errno_t get_rapidrate(double *rapid_rate);
352
360 errno_t set_tool_data(int id, const CartesianPose *tcp, const char *name);
361
367 errno_t set_tool_id(const int id);
368
374 errno_t get_tool_id(int *id);
375
382 errno_t get_tool_data(int id, CartesianPose *tcp);
383
391 errno_t set_user_frame_data(int id, const CartesianPose *user_frame, const char *name);
392
398 errno_t set_user_frame_id(const int id);
399
405 errno_t get_user_frame_id(int *id);
406
413 errno_t get_user_frame_data(int id, CartesianPose *tcp);
414
420 errno_t drag_mode_enable(BOOL enable);
421
427 errno_t is_in_drag_mode(BOOL *in_drag);
428
435
441 errno_t get_tcp_position(CartesianPose *tcp_position);
442
448 errno_t get_joint_position(JointValue *joint_position);
449
455 errno_t is_in_collision(BOOL *in_collision);
456
462 errno_t is_on_limit(BOOL *on_limit);
463
469 errno_t is_in_pos(BOOL *in_pos);
470
477 errno_t set_in_pos_thresholding(const double thresholding);
478
485 errno_t get_in_pos_thresholding(double *thresholding);
486
492
497 errno_t clear_error();
498
504 errno_t set_collision_level(const int level);
505
510 errno_t get_collision_level(int *level);
511
512 // /**
513 // * @brief
514 // * @param
515 // * @return ERR_SUCC 成功 其他失败
516 // */
517 // errno_t set_collision_option(CollisionOption option, CollisionOptionSettingType type = CollisionOptionSettingType::CollitionOption_ReboundAngle);
518
519
527 errno_t kine_inverse(const JointValue *ref_pos, const CartesianPose *cartesian_pose, JointValue *joint_pos);
528
535 errno_t kine_forward(const JointValue *joint_pos, CartesianPose *cartesian_pose);
536
543 errno_t rpy_to_rot_matrix(const Rpy *rpy, RotMatrix *rot_matrix);
544
551 errno_t rot_matrix_to_rpy(const RotMatrix *rot_matrix, Rpy *rpy);
552
559 errno_t quaternion_to_rot_matrix(const Quaternion *quaternion, RotMatrix *rot_matrix);
560
567 errno_t rot_matrix_to_quaternion(const RotMatrix *rot_matrix, Quaternion *quaternion);
568
574 errno_t set_error_handler(CallBackFuncType func);
575
581 errno_t set_payload(const PayLoad *payload);
582
588 errno_t get_payload(PayLoad *payload);
589
595 errno_t get_sdk_version(char *version);
596
603 errno_t get_controller_ip(char *controller_name, char *ip_list);
604
611
616 errno_t motion_abort();
617
622 errno_t set_errorcode_file_path(char *path);
623
628 errno_t get_last_error(ErrorCode *code);
629
634 errno_t set_debug_mode(BOOL mode);
635
641 errno_t set_traj_config(const TrajTrackPara *para);
642
649
656 errno_t set_traj_sample_mode(const BOOL mode, char *filename);
657
663 errno_t get_traj_sample_status(BOOL *sample_status);
664
671
678 errno_t rename_traj_file_name(const char *src, const char *dest);
679
685 errno_t remove_traj_file(const char *filename);
686
692 errno_t generate_traj_exe_file(const char *filename);
693
699
705 errno_t servo_move_use_joint_LPF(double cutoffFreq);
706
714 errno_t servo_move_use_joint_NLF(double max_vr, double max_ar, double max_jr);
715
726 errno_t servo_move_use_carte_NLF(double max_vp, double max_ap, double max_jp, double max_vr, double max_ar, double max_jr);
727
736 errno_t servo_move_use_joint_MMF(int max_buf, double kp, double kv, double ka);
737
744 errno_t servo_speed_foresight(int max_buf, double kp);
745
752 static errno_t static_Get_SDK_filepath(char* path, int size);
753
760 errno_t get_SDK_filepath(char* path, int size);
761
767 errno_t set_SDK_filepath(const char *filepath);
768
772 static errno_t static_Set_SDK_filepath(const char *filepath);
773
779 errno_t set_torsenosr_brand(int sensor_brand);
780
786 errno_t get_torsenosr_brand(int *sensor_brand);
787
793 errno_t set_torque_sensor_mode(int sensor_mode);
794
805 errno_t set_admit_ctrl_config(int axis, int opt, double ftUser, double ftConstant, int ftNnormalTrack, double ftReboundFK);
806
813
819 errno_t get_torq_sensor_identify_staus(int *identify_status);
820
827
833 errno_t set_torq_sensor_tool_payload(const PayLoad *payload);
834
841
847 errno_t enable_admittance_ctrl(const int enable_flag);
848
855 errno_t set_compliant_type(int sensor_compensation, int compliance_type);
856
863 errno_t get_compliant_type(int *sensor_compensation, int *compliance_type);
864
870 errno_t get_admit_ctrl_config(RobotAdmitCtrl *admit_ctrl_cfg);
871
879 errno_t set_torque_sensor_comm(const int type, const char *ip_addr, const int port);
880
888 errno_t get_torque_sensor_comm(int *type, char *ip_addr, int *port);
889
894 errno_t set_torque_sensor_filter(const float torque_sensor_filter);
895
900 errno_t get_torque_sensor_filter(float *torque_sensor_filter);
901
906 errno_t set_torque_sensor_soft_limit(const FTxyz torque_sensor_soft_limit);
907
912 errno_t get_torque_sensor_soft_limit(FTxyz *torque_sensor_soft_limit);
913
919
925 errno_t set_vel_compliant_ctrl(const VelCom *vel_cfg);
926
932 errno_t set_compliance_condition(const FTxyz *ft);
933
940 errno_t set_network_exception_handle(float millisecond, ProcessType mnt);
941
947 errno_t set_status_data_update_time_interval(float millisecond);
948
954 errno_t set_block_wait_timeout(float seconds);
955
961 errno_t set_ft_ctrl_frame(const int ftFrame);
962
968 errno_t get_ft_ctrl_frame(int* ftFrame);
969
975 errno_t get_dh_param(DHParam* dh_param);
976
983 errno_t set_installation_angle(double angleX, double angleZ);
984
991 errno_t get_installation_angle(Quaternion* quat, Rpy* appang);
992
999 errno_t set_tio_vout_param(int vout_enable, int vout_vol);
1000
1007 errno_t get_tio_vout_param(int* vout_enable, int* vout_vol);
1008
1014 errno_t add_tio_rs_signal(SignInfo sign_info);
1015
1021 errno_t del_tio_rs_signal(const char* sig_name);
1022
1029 errno_t send_tio_rs_command(int chn_id, uint8_t* data,int buffsize);
1030
1036 errno_t get_rs485_signal_info(SignInfo* sign_info_array, int* array_len);
1037
1046 errno_t set_tio_pin_mode(int pin_type, int pin_mode);
1047
1056 errno_t get_tio_pin_mode(int pin_type, int* pin_mode);
1057
1063 errno_t set_rs485_chn_comm(ModRtuComm mod_rtu_com);
1064
1070 errno_t get_rs485_chn_comm(ModRtuComm* mod_rtu_com);
1071
1078 errno_t set_rs485_chn_mode(int chn_id, int chn_mode);
1079
1086 errno_t get_rs485_chn_mode(int chn_id, int* chn_mode);
1087
1093
1099 errno_t init_ftp_client_with_ssl(char* password);
1100
1113 errno_t download_file(char* local, char* remote, int opt);
1114
1122 errno_t upload_file(char* local, char* remote, int opt);
1123
1124
1131 errno_t del_ftp_file(char* remote, int opt);
1132
1140 errno_t rename_ftp_file(char* remote, char* des, int opt);
1141
1149 errno_t get_ftp_dir(const char* remotedir, int type, char* ret);
1150
1151 ~JAKAZuRobot();
1152
1153
1154
1155private:
1156 class BIFClass;
1157 BIFClass *ptr;
1158};
1159
1160
1161#undef DLLEXPORT_API
1162#endif
Definition JAKAZuRobot.h:50
errno_t init_ftp_client_with_ssl(char *password)
与控制器建立加密ftp链接(需要app登录且控制器版本支持)
errno_t servo_p(const CartesianPose *cartesian_pose, MoveMode move_mode)
机器人笛卡尔空间位置控制模式
errno_t get_user_frame_data(int id, CartesianPose *tcp)
查询使用的用户坐标系信息
errno_t set_installation_angle(double angleX, double angleZ)
设置安装角度
errno_t get_ft_ctrl_frame(int *ftFrame)
获取导纳控制运动坐标系
errno_t get_loaded_program(char *file)
获取已加载的作业程序名字
errno_t power_off()
关闭机器人电源
errno_t login_out()
断开控制器连接
errno_t servo_speed_foresight(int max_buf, double kp)
SERVO模式下速度前瞻参数设置
errno_t get_installation_angle(Quaternion *quat, Rpy *appang)
获取安装角度
errno_t set_compliance_condition(const FTxyz *ft)
设置柔顺控制力矩条件
errno_t get_last_error(ErrorCode *code)
获取机器人运行过程中最后一个错误码,当调用clear_error时,最后一个错误码会清零
errno_t get_program_state(ProgramState *status)
获取机器人作业程序执行状态
errno_t disable_force_control()
关闭力控
errno_t program_pause()
暂停当前运行的作业程序
errno_t program_abort()
终止当前执行的作业程序
errno_t servo_move_use_none_filter()
SERVO模式下不使用滤波器,该指令在SERVO模式下不可设置,退出SERVO后可设置
errno_t shut_down()
机器人控制柜关机
errno_t servo_j(const JointValue *joint_pos, MoveMode move_mode)
机器人关节空间位置控制模式
errno_t get_sdk_version(char *version)
获取SDK版本号
errno_t rpy_to_rot_matrix(const Rpy *rpy, RotMatrix *rot_matrix)
欧拉角到旋转矩阵的转换
errno_t rot_matrix_to_rpy(const RotMatrix *rot_matrix, Rpy *rpy)
旋转矩阵到欧拉角的转换
errno_t set_digital_output(IOType type, int index, BOOL value)
设置数字输出变量(DO)的值
errno_t get_current_line(int *curr_line)
获取当前机器人作业程序的执行行号
errno_t rename_traj_file_name(const char *src, const char *dest)
重命名轨迹复现数据的文件名
errno_t set_rapidrate(double rapid_rate)
设置机器人运行倍率
errno_t get_torque_sensor_soft_limit(FTxyz *torque_sensor_soft_limit)
获取力传感器的传感器限位参数配置
errno_t disable_robot()
控制机器人下使能
errno_t servo_move_use_joint_NLF(double max_vr, double max_ar, double max_jr)
SERVO模式下关节空间非线性滤波,该指令在SERVO模式下不可设置,退出SERVO后可设置
errno_t set_torque_sensor_mode(int sensor_mode)
开启或关闭力矩传感器
errno_t set_ft_ctrl_frame(const int ftFrame)
设置导纳控制运动坐标系
errno_t set_payload(const PayLoad *payload)
机器人负载设置
errno_t set_in_pos_thresholding(const double thresholding)
设置机器人运动判断inpos的阈值,默认为0.003rad
errno_t set_user_frame_id(const int id)
设置当前使用的用户坐标系ID
errno_t close_ftp_client()
断开与控制器ftp链接
errno_t servo_p(const CartesianPose *cartesian_pose, MoveMode move_mode, unsigned int step_num)
机器人笛卡尔空间位置控制模式
errno_t kine_forward(const JointValue *joint_pos, CartesianPose *cartesian_pose)
计算指定关节位置在当前工具、当前安装角度以及当前用户坐标系设置下的位姿值
errno_t get_tool_data(int id, CartesianPose *tcp)
查询使用的工具信息
errno_t upload_file(char *local, char *remote, int opt)
从控制器上传指定类型和名称的文件到本地
errno_t servo_move_use_joint_MMF(int max_buf, double kp, double kv, double ka)
SERVO模式下关节空间多阶均值滤波器,该指令在SERVO模式下不可设置,退出SERVO后可设置
errno_t get_torque_sensor_comm(int *type, char *ip_addr, int *port)
获取力控传感器ip地址
errno_t kine_inverse(const JointValue *ref_pos, const CartesianPose *cartesian_pose, JointValue *joint_pos)
计算指定位姿在当前工具、当前安装角度以及当前用户坐标系设置下的逆解
errno_t get_rs485_chn_comm(ModRtuComm *mod_rtu_com)
RS485通讯参数查询
errno_t get_tio_pin_mode(int pin_type, int *pin_mode)
获取tio模式
errno_t set_torsenosr_brand(int sensor_brand)
设置传感器品牌
errno_t get_tcp_position(CartesianPose *tcp_position)
获取当前设置下工具末端的位姿
errno_t program_resume()
继续运行当前暂停的作业程序
errno_t program_run()
运行当前加载的作业程序
errno_t servo_move_use_carte_NLF(double max_vp, double max_ap, double max_jp, double max_vr, double max_ar, double max_jr)
SERVO模式下笛卡尔空间非线性滤波,该指令在SERVO模式下不可设置,退出SERVO后可设置
errno_t get_compliant_type(int *sensor_compensation, int *compliance_type)
获取力控类型和传感器初始化状态
errno_t set_user_frame_data(int id, const CartesianPose *user_frame, const char *name)
设置指定编号的用户坐标系信息
errno_t get_joint_position(JointValue *joint_position)
获取当前机器人关节角度
errno_t generate_traj_exe_file(const char *filename)
控制器中轨迹复现数据文件生成控制器执行脚本
errno_t get_exist_traj_file_name(MultStrStorType *filename)
查询控制器中已经存在的轨迹复现数据的文件名
errno_t set_torq_sensor_tool_payload(const PayLoad *payload)
设置传感器末端负载
errno_t is_extio_running(BOOL *is_running)
查询扩展IO模块是否运行
errno_t get_SDK_filepath(char *path, int size)
get SDK log path
errno_t set_torque_sensor_filter(const float torque_sensor_filter)
设置力控的低通滤波器的值
errno_t joint_move(const JointValue *joint_pos, MoveMode move_mode, BOOL is_block, double speed)
机器人关节运动
errno_t set_tio_vout_param(int vout_enable, int vout_vol)
设置tioV3电压参数
errno_t set_tool_id(const int id)
设置当前使用的工具ID
errno_t remove_traj_file(const char *filename)
删除控制器中轨迹复现数据文件
errno_t get_controller_ip(char *controller_name, char *ip_list)
获取控制器IP
errno_t rot_matrix_to_quaternion(const RotMatrix *rot_matrix, Quaternion *quaternion)
旋转矩阵到四元数的转换
errno_t get_rapidrate(double *rapid_rate)
获取机器人运行倍率
errno_t set_errorcode_file_path(char *path)
设置错误码文件路径,需要使用get_last_error接口时需要设置错误码文件路径,如果不使用get_last_error接口,则不需要设置该接口
errno_t get_rs485_chn_mode(int chn_id, int *chn_mode)
RS485通讯模式查询
errno_t start_torq_sensor_payload_identify(const JointValue *joint_pos)
开始辨识工具末端负载
errno_t get_tio_vout_param(int *vout_enable, int *vout_vol)
获取tioV3电压参数
errno_t get_analog_input(IOType type, int index, float *result)
获取模拟量输入变量(AI)的值
errno_t init_ftp_client()
与控制器建立ftp链接
errno_t add_tio_rs_signal(SignInfo sign_info)
添加或修改信号量
errno_t set_admit_ctrl_config(int axis, int opt, double ftUser, double ftConstant, int ftNnormalTrack, double ftReboundFK)
设置柔顺控制参数
errno_t get_analog_output(IOType type, int index, float *result)
获取模拟量输出变量(AO)的值
errno_t set_traj_sample_mode(const BOOL mode, char *filename)
采集轨迹复现数据控制开关
static errno_t static_Get_SDK_filepath(char *path, int size)
get SDK log path
errno_t clear_error()
错误状态清除
errno_t is_in_drag_mode(BOOL *in_drag)
查询机器人是否处于拖拽模式
errno_t rename_ftp_file(char *remote, char *des, int opt)
重命名控制器指定类型和名称的文件
errno_t linear_move(const CartesianPose *end_pos, MoveMode move_mode, BOOL is_block, double speed, double accel, double tol, const OptionalCond *option_cond, double ori_vel=3.14, double ori_acc=12.56)
机器人末端直线运动
errno_t get_rs485_signal_info(SignInfo *sign_info_array, int *array_len)
获取信号量信息
errno_t get_traj_config(TrajTrackPara *para)
获取轨迹复现配置参数
errno_t program_load(const char *file)
加载指定的作业程序
errno_t del_tio_rs_signal(const char *sig_name)
删除信号量
errno_t get_user_frame_id(int *id)
查询当前使用的用户坐标系ID
errno_t set_status_data_update_time_interval(float millisecond)
设置机器人状态数据自动更新时间间隔
errno_t get_traj_sample_status(BOOL *sample_status)
采集轨迹复现数据状态查询
errno_t get_robot_state(RobotState *state)
获取机器人状态
errno_t get_admit_ctrl_config(RobotAdmitCtrl *admit_ctrl_cfg)
获取力控柔顺控制参数
errno_t jog(int aj_num, MoveMode move_mode, CoordType coord_type, double vel_cmd, double pos_cmd)
控制机器人手动模式下运动
errno_t drag_mode_enable(BOOL enable)
控制机器人进入或退出拖拽模式
errno_t servo_j(const JointValue *joint_pos, MoveMode move_mode, unsigned int step_num)
机器人关节空间位置控制模式
errno_t enable_admittance_ctrl(const int enable_flag)
力控拖拽使能
errno_t get_digital_input(IOType type, int index, BOOL *result)
查询数字输入(DI)状态
errno_t get_robot_status(RobotStatus *status)
获取机器人状态数据
errno_t set_network_exception_handle(float millisecond, ProcessType mnt)
设置网络异常,SDK与机器人控制器失去连接后多长时间机器人控制器终止机械臂当前运动
errno_t get_tool_id(int *id)
查询当前使用的工具ID
errno_t quaternion_to_rot_matrix(const Quaternion *quaternion, RotMatrix *rot_matrix)
四元数到旋转矩阵的转换
errno_t collision_recover()
碰撞之后从碰撞保护模式恢复
errno_t get_dh_param(DHParam *dh_param)
获取dh参数
errno_t set_error_handler(CallBackFuncType func)
注册机器人出现错误时的回调函数
errno_t set_tio_pin_mode(int pin_type, int pin_mode)
设置tio模式
errno_t servo_move_use_joint_LPF(double cutoffFreq)
SERVO模式下关节空间一阶低通滤波,该指令在SERVO模式下不可设置,退出SERVO后可设置
errno_t set_debug_mode(BOOL mode)
设置是否开启调试模式,选择TRUE时,开始调试模式,此时会在标准输出流中输出调试信息,选择FALSE时,不输出调试信息
errno_t set_torque_sensor_comm(const int type, const char *ip_addr, const int port)
设置力控传感器ip地址
errno_t power_on()
errno_t servo_move_enable(BOOL enable)
机器人SERVO MOVE模式使能
errno_t get_collision_level(int *level)
获取机器人设置的碰撞等级
errno_t set_traj_config(const TrajTrackPara *para)
设置轨迹复现配置参数
errno_t joint_move(const JointValue *joint_pos, MoveMode move_mode, BOOL is_block, double speed, double acc, double tol, const OptionalCond *option_cond)
机器人关节运动
errno_t del_ftp_file(char *remote, int opt)
从控制器删除指定类型和名称的文件
errno_t get_in_pos_thresholding(double *thresholding)
获取机器人运动判断inpos的阈值,默认为0.003rad
errno_t linear_move(const CartesianPose *end_pos, MoveMode move_mode, BOOL is_block, double speed)
机器人末端直线运动
errno_t is_in_pos(BOOL *in_pos)
查询机器人运动是否停止
errno_t login_in(const char *ip)
创建机器人控制句柄
errno_t set_collision_level(const int level)
设置机器人碰撞等级
errno_t motion_abort()
终止当前机械臂运动
errno_t get_torq_sensor_payload_identify_result(PayLoad *payload)
获取末端负载辨识结果
errno_t set_rs485_chn_mode(int chn_id, int chn_mode)
RS485通讯模式配置
errno_t send_tio_rs_command(int chn_id, uint8_t *data, int buffsize)
RS485发送命令
errno_t get_torsenosr_brand(int *sensor_brand)
获取传感器品牌
errno_t jog_stop(int num)
控制机器人手动模式下运动停止
errno_t set_torque_sensor_soft_limit(const FTxyz torque_sensor_soft_limit)
设置力传感器的传感器限位参数配置
errno_t get_torq_sensor_tool_payload(PayLoad *payload)
获取传感器末端负载
errno_t set_vel_compliant_ctrl(const VelCom *vel_cfg)
设置速度柔顺控制参数
errno_t set_analog_output(IOType type, int index, float value)
设置模拟输出变量的值(AO)的值
JAKAZuRobot()
机械臂控制类构造函数
errno_t get_torq_sensor_identify_staus(int *identify_status)
获取末端负载辨识状态
errno_t set_tool_data(int id, const CartesianPose *tcp, const char *name)
设置指定编号的工具信息
errno_t circular_move(const CartesianPose *end_pos, const CartesianPose *mid_pos, MoveMode move_mode, BOOL is_block, double speed, double accel, double tol, const OptionalCond *option_cond, int circle_cnt=0, int circle_mode=0)
机器人末端圆弧运动
errno_t get_torque_sensor_filter(float *torque_sensor_filter)
获取力控的低通滤波器的值
errno_t download_file(char *local, char *remote, int opt)
从控制器下载指定类型和名称的文件到本地
errno_t get_digital_output(IOType type, int index, BOOL *result)
查询数字输出(DO)状态
errno_t is_on_limit(BOOL *on_limit)
查询机器人是否超出限位
errno_t get_ftp_dir(const char *remotedir, int type, char *ret)
查询控制器目录
errno_t enable_robot()
控制机器人上使能
errno_t is_in_collision(BOOL *in_collision)
查询机器人是否处于碰撞保护模式
errno_t set_rs485_chn_comm(ModRtuComm mod_rtu_com)
RS485通讯参数配置
errno_t set_block_wait_timeout(float seconds)
设置机器人阻塞等待超时时间
static errno_t static_Set_SDK_filepath(const char *filepath)
同set_SDK_filepath
errno_t set_SDK_filepath(const char *filepath)
设置SDK日志路径
errno_t set_compliant_type(int sensor_compensation, int compliance_type)
设置力控类型和传感器初始化状态
errno_t get_payload(PayLoad *payload)
获取机器人负载数据
笛卡尔空间位姿类型
Definition jktypes.h:52
DH参数
Definition jktypes.h:377
机器人错误码数据类型
Definition jktypes.h:271
力传感器的受力分量和力矩分量
Definition jktypes.h:355
关节位置数据类型
Definition jktypes.h:125
rs485RTU配置参数
Definition jktypes.h:401
多个字符串存储数据类型
Definition jktypes.h:292
运动参数可选项
Definition jktypes.h:301
负载数据类型
Definition jktypes.h:116
四元数姿态数据类型
Definition jktypes.h:41
机器人柔顺控制参数类型
Definition jktypes.h:331
机器人状态数据
Definition jktypes.h:166
机器人状态监测数据,使用get_robot_status函数更新机器人状态数据
Definition jktypes.h:236
旋转矩阵数据类型
Definition jktypes.h:61
欧拉角姿态数据类型
Definition jktypes.h:31
rs485信号量参数
Definition jktypes.h:388
轨迹复现配置参数存储数据类型
Definition jktypes.h:280
速度柔顺控制等级和比率等级设置 速度柔顺控制分三个等级,并且 1>rate1>rate2>rate3>rate4>0 等级为1时,只能设置rate1,rate2两个等级。rate3,...
Definition jktypes.h:343